Skip to content


ai  101  pytorch  classification  nvidia  cuda  install  tensorrt  yolo  ardupilot  None  ros2  dds  micro ros  xrce  sitl  plugin  SITL  debug  rangefinder  pymavlink  mavros  gazebo  distance sensor  system_time  timesync  cmake  gtest  ctest  cpp  c++  format  fmt  multithreading  spdlog  camera  coordinate system  orb  matching  opencv  build  transformation  computer vision  homography  optical flow  of  trackers  cv  cyclonedds  eprosima  fastdds  simulation  config  ignition  bridge  sdf  tips  ign-transport  sensors  lidar  aptly  apt  encryption  pgp  docker  git  bundle  github  hooks  pre-commit  lxd  container  lxc  x11  profile  vscode  marpit  presentation  marp  markdown  mermaid  video  ffmpeg  gstreamer  cheat-sheet  sdp  v4l2loopback  gi  snippets  cheat Sheet  python  asyncio  future  click  cli  numpy  project  template  black  isort  docs  project document  docstrings  flake8  linter  git-hook  mypy  unittest  pytest  pylint  mock  iterator  generator  logging  tuple  namedtuple  typing  annotation  pyzmq  zmq  msgpack  action  namespace  remap  control2  ros2_control  gdb  qos  tag  plugins  msg  node  zero-copy  shm  tutorial  algorithm  calibration  diff  pid  dev  colcon  colcon_cd  rpi  arm  qemu  settings  behavior  plot  visualization  debugging  diagnostic  diagnostics  tutorials  gst  math  apm  rat_runtime_monitor  web  rosbridge  vue  binding  discovery  gazebo-classic  launch  spawn  cook  gps  imu  ray  gazebo_ros_ray_sensor  ultrsonic  range  ultrasonic  gazebo classic  wrench  effort  odom  ign  gz  xacro  ros_ign  diff_drive  odometry  joint_state  argument  OpaqueFunction  DeclareLaunchArgument  LaunchConfiguration  tmux  nav  slam  test  rclpy  executor  MultiThreadedExecutor  SingleThreadedExecutor  param  dynamic-reconfigure  service  client  setup.py  package.xml  parameter  parameters  custom  msgs  executers  pub  sub  rqt  rviz  rviz2  pose  marker  tf2  deb  package  setup  local_setup  rosdep  package manager  project settings  vcstool  cross-compiler  nano  texture  tmuxp  rootfs  embedded  zah  linux  rm  ubuntu  ip  ss  network  netstat  snap  deploy  ssh  systemd  mkdocs  extensions  socat  networking  serial  udp  tc  mtu  select  px4  robotics  kalman_filter  kalman  filter  control  todo  vscode-ext  json  yaml  schema  yocto  poky  world  gazebo_ros2_control  position_controller  effort_controller  velocity_controller  urdf  gazebo_ros_force  gazebo_ros_joint_state_publisher  robot_state_publisher  joint_state_publisher  projects  vrx  buoyancy 

ROS2 Params node control


ParameterDescriptor#

Code#

  • Add parameter descriptor
    • Add range validator
  • Add add_on_set_parameter_callback
param_control.py
import rclpy
from rclpy.node import Node
from rcl_interfaces.msg import SetParametersResult
from rcl_interfaces.msg import ParameterDescriptor, IntegerRange, ParameterType
from rclpy.parameter import Parameter
from typing import List

class BasicParams(Node):
    def __init__(self):
        super().__init__('basic_param')
        self.get_logger().info("param control")

        my_int_descriptor = ParameterDescriptor(
            description="my int param",
            type=ParameterType.PARAMETER_INTEGER
        )
        range = IntegerRange(from_value=10, to_value=110)
        my_int_descriptor.integer_range.append(range)
        self.declare_parameter('my_int', value=100, descriptor=my_int_descriptor)

        self.my_int = self.get_parameter("my_int").value

        self.add_on_set_parameters_callback(self.__parameters_handler)

    def __parameters_handler(self, params: List[Parameter]):
        success = True
        for param in params:
            self.get_logger().info(param.name)
            self.get_logger().info(str(param.value))
        return SetParametersResult(successful=success)

def main(args=None):
    rclpy.init(args=args)
    node = BasicParams()
    rclpy.spin(node)
    node.destroy_node()
    rclpy.shutdown()

if __name__ == "__main__":
    main()

usage#

ros2 param set /basic_param my_int 100
#
Set parameter successful

ros2 param set /basic_param my_int 120
#
Setting parameter failed: Parameter my_int out of range. Min: 10, Max: 110, value: 120

ros2 param set /basic_param my_int 1
#
Setting parameter failed: Parameter my_int out of range. Min: 10, Max: 110, value: 1

rqt_reconfigure#

ros2 run rqt_reconfigure rqt_reconfigure


add_on_set_parameters_callback#

The function that is called whenever parameters are set for the node

Demo#

Using add_on_set_parameters_callback to run validation

import rclpy
from rclpy.node import Node
from rcl_interfaces.msg import SetParametersResult
from rcl_interfaces.msg import ParameterDescriptor, IntegerRange, ParameterType
from rclpy.parameter import Parameter
from typing import List

class BasicParams(Node):
    def __init__(self):
        super().__init__('basic_param')
        self.get_logger().info("param control")

        my_int_descriptor = ParameterDescriptor(
            description="my int param",
            type=ParameterType.PARAMETER_INTEGER
        )

        self.declare_parameter('my_int', value=100, descriptor=my_int_descriptor)

        self.my_int = self.get_parameter("my_int").value


        self.add_on_set_parameters_callback(self.__parameters_handler)

    def __parameters_handler(self, params: List[Parameter]):
        success = True
        for param in params:
            if param.name == "my_int":
                if param.value > 50:
                    success = False
        return SetParametersResult(successful=success)

def main(args=None):
    rclpy.init(args=args)
    node = BasicParams()
    rclpy.spin(node)
    node.destroy_node()
    rclpy.shutdown()

if __name__ == "__main__":
    main()

usage#

# Set successful
ros2 param set /basic_param my_int 1
Set parameter successful

# Set Failed
ros2 param set /basic_param my_int 100
Setting parameter failed

# Read again
ros2 param get /basic_param my_int
Integer value is: 1

rqt_reconfigure#

ros2 run rqt_reconfigure rqt_reconfigure